Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix map display for moving TF frame #483

Merged
merged 1 commit into from
Dec 2, 2019
Merged

Fix map display for moving TF frame #483

merged 1 commit into from
Dec 2, 2019

Conversation

jacobperron
Copy link
Member

Instead of the current time, use Time(0) to get the latest available transform as a fallback.
This is the same logic that is applied in RViz from ROS 1.

Resolves #332

Although we are using TF message_filters to deliver the map to the display, the display itself is doing a transformation:

if (!context_->getFrameManager()->transform(frame_, transform_time, current_map_.info.origin,
position, orientation) &&
!context_->getFrameManager()->transform(frame_, context_->getClock()->now(),
current_map_.info.origin, position, orientation))

And even though it is using the current time (just a few lines before), it is off by less than a second causing the extrapolation exception. I noticed the ROS 1 implementation is slightly different, defaulting to the latest available transform by passing Time(0) (the related PR is ros-visualization/rviz#1066):

  if (!context_->getFrameManager()->transform(frame_, transform_time, current_map_.info.origin, position, orientation) &&
      !context_->getFrameManager()->transform(frame_, ros::Time(0), current_map_.info.origin, position, orientation))

https://github.com/ayrton04/rviz/blob/8f482f494ee4031ed04b3065a9755710b61176bf/src/rviz/default_plugin/map_display.cpp#L719-L720

Instead of the current time, use Time(0) to get the latest available transform as a fallback.
This is the same logic that is applied in RViz from ROS 1.

Resolves #332

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
@jacobperron
Copy link
Member Author

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

@jacobperron
Copy link
Member Author

IT'S ALIVE!
rviz_332

@jacobperron jacobperron added the in review Waiting for review (Kanban column) label Nov 27, 2019
@Martin-Idel
Copy link
Contributor

I guess using Time(0) should be the same in all displays? If that is true, a quick search reveals that this is also wrong in the axes display (my bad) and all pointcloud displays (see pointcloud common). The background is that when we ported most of the displays, the time API wasn't finished and we mostly tested with static publishers.

Should this be done in a different ticket or do you prefer to do it here?

@jacobperron
Copy link
Member Author

Should this be done in a different ticket or do you prefer to do it here?

I also noticed these other occurrences. I was going to investigate further to see if I can reproduce the same issue with the other displays before proceeding. I can create a ticket for (potentially) fixing the other displays.

@jacobperron
Copy link
Member Author

I've opened up a follow-up #484

Copy link
Member

@wjwwood wjwwood left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

lgtm, thanks for looking into it!

@wjwwood wjwwood merged commit d95bf16 into ros2 Dec 2, 2019
@wjwwood wjwwood deleted the jacob/fix_332 branch December 2, 2019 20:56
jacobperron added a commit that referenced this pull request Jul 20, 2020
Instead of the current time, use Time(0) to get the latest available transform as a fallback.
This is the same logic that is applied in RViz from ROS 1.

Resolves #332

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
jacobperron added a commit that referenced this pull request Jul 20, 2020
Instead of the current time, use Time(0) to get the latest available transform as a fallback.
This is the same logic that is applied in RViz from ROS 1.

Resolves #332

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
jacobperron added a commit that referenced this pull request Jul 22, 2020
Instead of the current time, use Time(0) to get the latest available transform as a fallback.
This is the same logic that is applied in RViz from ROS 1.

Resolves #332

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
jacobperron added a commit that referenced this pull request Oct 27, 2020
Instead of the current time, use Time(0) to get the latest available transform as a fallback.
This is the same logic that is applied in RViz from ROS 1.

Resolves #332

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
in review Waiting for review (Kanban column)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

laser scans not showing when fixed frame is not equal to the laser scans frame id
3 participants